(!) Please ask about problems and questions regarding this tutorial on answers.ros.org. Don't forget to include in your question the link to this page, the versions of your OS & ROS, and also add appropriate tags.

Loading and detecting previously learned templates

Description: In this tutorial we learn how to write a program that loads and detects templates.

Tutorial Level: BEGINNER

Overall structure

For this task we use three nodes, the one which we will write in the following (and which is already available in fast_template_detector/src/detectors/multi_class_candidate_detector.cpp), the gradient_discretizer (see fast_template_detector/src/discretizers/gradient_discretizer.cpp) and the candidate_visualizer (see fast_template_detector/src/visualizers/candidate_visualizer.cpp).

The gradient_discretizer

The gradient_discretizer subscribes for an image (/narrow_stereo/left/image_raw by default if the script fast_template_detector/run_gradient_discretize.sh is used to run it) and publishes a DiscretizedData message for each image which contains the binary data.

The detector

The detector will subscribe for DiscretizedData, which is used for detecting the learned templates. The detected instances of the stored templates are published in a DetectionCandidates message.

The candidate_visualizer

The candidate_visualizer subscribes for an image and for DetectionCandidates. The detected instances supplied by the DetectionCandidates message are simply visualized in the corresponding image.

The code

In the following we explain the code of the learner which can be found in fast_template_detector/src/detectors/multi_class_candidate_detector.cpp. In the following we discuss the single parts of it.

The main function

int
main(
  int argc,
  char ** argv )
{
  cvNamedWindow ( "Image Window", CV_WINDOW_AUTOSIZE );

  ::ros::init (argc, argv, "multi_class_candidate_detector");
  ::ros::NodeHandle nodeHandle;
  
  MultiClassCandidateDetector detector (
    nodeHandle, 
    (argc > 1) ? argv[1] : "test.ftd", 
    (argc > 2) ? atoi (argv[2]) : 80, 
    (argc > 3) ? argv[3] : "raw");
  
  ::ros::spin ();
}

In the main function we first initialize the ros system and create a new node handle. Then we create the detector, where we specify the name of the file used to load the stored templates and the threshold used to decide whether a template is detected at a certain position. The threshold specifies the percentage (0-100) of the maximum possible matching response.

The constructor

class MultiClassCandidateDetector
{

public:
  
  MultiClassCandidateDetector (
    ros::NodeHandle & nh,
    const std::string& templateFileName, 
    const int threshold,
    const std::string& transport )
  {
    std::string topic = nh.resolveName("discretized_data");
  
    dataSubscriber_ = nh.subscribe<fast_template_detector::DiscretizedData> (
      topic, 1, &MultiClassCandidateDetector::detect, this);
    candidatePublisher_ = nh.advertise<fast_template_detector::DetectionCandidates> (
      "detection_candidates", 100);
    
    threshold_ = threshold;
    
    const int regionSize = 7;
    const int templateHorizontalSamples = 154/regionSize;
    const int templateVerticalSamples = 154/regionSize;
    const int numOfCharsPerElement = 1;
    
    templateDetector_ = new ::ftd::FastTemplateDetectorVS (
      templateHorizontalSamples, 
      templateVerticalSamples, 
      regionSize, 
      numOfCharsPerElement, 
      10);
    
    templateDetector_->load(templateFileName);
  }
  
  ~MultiClassCandidateDetector ()
  {
    delete templateDetector_;
  }

private:

  int threshold_;

  ::ros::Subscriber dataSubscriber_;
  ::ros::Publisher candidatePublisher_;
  ::sensor_msgs::CvBridge bridge_;
  
  ::ftd::FastTemplateDetectorVS * templateDetector_;
  
};

In the constructor we first setup the subscriber for the DiscretizedData and the publisher for the DetectionCandidates. Then we specify the size of the template and the size of each discretization bin and use this information to setup the template detector. After this, we load the stored templates.

The detect function

  void 
    detect(
      const ::fast_template_detector::DiscretizedDataConstPtr & dataMsg )
  {
    ROS_INFO("Received data"); 
        
    // copy data
    const int horizontalSamples = dataMsg->horizontalSamples;
    const int verticalSamples = dataMsg->verticalSamples;
    const int regionWidth = dataMsg->binWidth;
    const int regionHeight = dataMsg->binHeight;
    
    unsigned char * data = new unsigned char[horizontalSamples*verticalSamples];
    
    int elementIndex = 0;
    for (std::vector<unsigned char>::const_iterator iter = dataMsg->data.begin (); 
    iter != dataMsg->data.end (); 
    ++iter)
    {
      data[elementIndex] = *iter;
      
      ++elementIndex;
    }
    
    // detect templates
    const int threshold = threshold_;
    
    const bool detectOnlyBestCandidatesPerPosition = false;
    std::list< ::ftd::Candidate* > * candidateList = templateDetector_->process(data, threshold, dataMsg->horizontalSamples, dataMsg->verticalSamples, detectOnlyBestCandidatesPerPosition);

    ::fast_template_detector::DetectionCandidates detectionCandidates;
    detectionCandidates.header.stamp = dataMsg->header.stamp;

    if (candidateList != NULL)
    {    
      for (int classIndex = 0; classIndex < templateDetector_->getNumOfClasses(); ++classIndex)
      {                 
        for (std::list< ::ftd::Candidate* >::iterator candidateIter = candidateList[classIndex].begin(); 
          candidateIter != candidateList[classIndex].end(); 
          ++candidateIter)
        {
          const int regionStartX = (*candidateIter)->getCol ();
          const int regionStartY = (*candidateIter)->getRow ();
                                                      
          ::fast_template_detector::DetectionCandidate candidate;
          candidate.response = (*candidateIter)->getMatchingResponse ();
          candidate.classId = classIndex;
          candidate.templateId = (*candidateIter)->getIndex ()-1;
          candidate.center.x = regionStartX+templateDetector_->getTemplateWidth ()/2;
          candidate.center.y = regionStartY+templateDetector_->getTemplateHeight ()/2;
          candidate.width = templateDetector_->getTemplateWidth ();
          candidate.height = templateDetector_->getTemplateHeight ();
            
          detectionCandidates.candidates.push_back (candidate);
        }
      }
                        
      for (int classIndex = 0; 
        classIndex < templateDetector_->getNumOfClasses(); 
        ++classIndex)
      {
        ::ftd::emptyPointerList(candidateList[classIndex]);
      }
      
      delete[] candidateList;
    }

    candidatePublisher_.publish(detectionCandidates);
    
    delete[] data;
  }

In the detect function we first copy the received data into an unsigned char array and pass this then to the detector. From this the detector returns a list of detection candidates. From these candidates we create the DetectionCandidates message to publish.

Compiling and Running the program

As stated before the source code of the presented program is already available in the SVN (see fast_template_detector/src/detectors/multi_class_candidate_detector.cpp). Therefore you only have to go to the fast_template_detector directory and run 'rosmake' to compile it:

$ rosmake

To run the program we need three consoles. In the first one we have to run the discretizer, e.g. a gradient discretizer:

$ ./run_gradient_discretizer.sh

In the second console we run the detector:

$ ./run_multi_class_candidate_detector.sh

And in the third one we run the visualizer:

$ ./run_candidate_visualizer.sh

The above scripts use the image data published as '/narrow_stereo/left/image_raw' for processing. If you want to use different image data you have to change the scripts.

Wiki: fast_template_detector/Tutorials/Loading and detecting previously saved templates (last edited 2010-08-24 08:21:31 by StefanHolzer)